9、RTAB-Map 3D mapping navigation

wiki:http://wiki.ros.org/rtabmap_ros

9.1、Introduction

This software package is the ROS function package of RTAB Map, which is an RGB-D SLAM method based on a global loop closure detector with real-time constraints. The software package can be used to generate a three-dimensional point cloud of the environment and create a two-dimensional occupancy grid map for navigation.

Overview

 

Start the command of the bottom layer, map building or navigation

lidar_type parameter: the type of lidar used: [a1, a2, a3, s1, s2].

Note: Astra + laser + Transbot is the fusion of depth camera and lidar; Astra + Transbot refers to pure vision, mainly using the function package depthimage_to_laserscan to convert the depth image into lidar data (the scanning range is different from lidar), and its mapping function Same as lidar.

Start visualization

View tf tree

Viewn node

Keyboard control node

9.2、Navigation

After starting up according to the above method, you can choose any method to control the map creation (handle control is recommended); the slower the map creation, the better the effect (especially the angular speed); the robot is full of the area to be created.

image-20210927112404927

When the map is completed, directly ctrl+c to exit the map node, the system will automatically save the map.

The default save path of the map is [~/.ros/rtabmap.db].

9.3、Navigation obstacle avoidance

Note: [R2] on the handle can cancel the target point.

When the navigation mode is turned on, the system automatically loads a 2D raster map, and cannot directly load a 3D map. It needs to be loaded manually.

image-20210927115122827

Load the 3D map (1, 2, 3), 4 is to add the rviz debugging tool.

image-20210927115230838

Steps for usage

9.4、Node rtabmap

9.4.1、Subscribed Topics

NameTypeAnalyze
odomnav_msgs/OdometryOdometry stream. Required if parameters subscribe_depth or subscribe_stereo are true and odom_frame_id is not set.
rgb/imagesensor_msgs/ImageRGB/Mono image
rgb/camera_infosensor_msgs/CameraInfoRGB camera metadata.
depth/imagesensor_msgs/ImageRegistered depth image.
scansensor_msgs/LaserScanLaser scan stream.
scan_cloudsensor_msgs/PointCloud2Laser scan point cloud stream.
left/image_rectsensor_msgs/ImageLeft RGB/Mono rectified image.
left/camera_infosensor_msgs/CameraInfoLeft camera metadata
right/image_rectsensor_msgs/ImageRight Mono rectified image.
right/camera_infosensor_msgs/CameraInfoRight camera metadata
goalgeometry_msgs/PoseStampedPlan a path to reach this goal using the current online map.
rgbd_imagertabmap_ros/RGBDImageRGB-D synchronized image, only when subscribe_rgbd is true.

9.4.2、Published Topics

NameTypeAnalyze
infortabmap_ros/InfoRTAB-Map's info.
mapDatartabmap_ros/MapDataRTAB-Map's graph and latest node data.
mapGraphrtabmap_ros/MapGraphRTAB-Map's graph only.
grid_mapnav_msgs/OccupancyGridOccupancy grid generated with laser scans
proj_mapnav_msgs/OccupancyGridDEPRECATED: use /grid_map topic instead with Grid/FromDepth=true.
cloud_mapsensor_msgs/PointCloud23D point cloud generated from the assembled local grids
cloud_obstaclessensor_msgs/PointCloud23D point cloud of obstacles generated from the assembled local grids
cloud_groundsensor_msgs/PointCloud23D point cloud of ground generated from the assembled local grids.
scan_mapsensor_msgs/PointCloud23D point cloud generated with the 2D scans or 3D scans
labelsvisualization_msgs/MarkerArrayConvenient way to show graph's labels in RVIZ.
global_pathnav_msgs/PathPoses of the planned global path. Published only once for each path planned.
local_pathnav_msgs/PathUpcoming local poses corresponding to those of the global path. Published on every map update.
goal_reachedstd_msgs/BoolStatus message if the goal is successfully reached or not.
goal_outgeometry_msgs/PoseStampedCurrent metric goal sent from the rtabmap's topological planner. For example, this can be connected move_base_simple/goal to move_base。
octomap_fulloctomap_msgs/OctomapGet an OctoMap. Available only if rtabmap_ros is built with octomap.
octomap_binaryoctomap_msgs/OctomapGet an OctoMap. Available only if rtabmap_ros is built with octomap.
octomap_occupied_spacesensor_msgs/PointCloud2A point cloud of the occupied space (obstacles and ground) of the OctoMap. Available only if rtabmap_ros is built with octomap.
octomap_obstaclessensor_msgs/PointCloud2A point cloud of the obstacles of the OctoMap. Available only if rtabmap_ros is built with octomap.
octomap_groundsensor_msgs/PointCloud2A point cloud of the ground of the OctoMap. Available only if rtabmap_ros is built with octomap.
octomap_empty_spacesensor_msgs/PointCloud2A point cloud of empty space of the OctoMap. Available only if rtabmap_ros is built with octomap.
octomap_gridnav_msgs/OccupancyGridThe projection of the OctoMap into a 2D occupancy grid map. Available only if rtabmap_ros is built with octomap.

9.4.3、Services

NameTypeAnalyze
get_maprtabmap_ros/GetMapCall this service to get the standard 2D occupancy grid
get_map_datartabmap_ros/GetMapCall this service to get the map data
publish_maprtabmap_ros/PublishMapCall this service to publish the map data
list_labelsrtabmap_ros/ListLabelsGet current labels of the graph.
update_parametersstd_srvs/EmptyThe node will update with current parameters of the rosparam server
resetstd_srvs/EmptyDelete the map
pausestd_srvs/EmptyPause mapping
resumestd_srvs/EmptyResume mapping
trigger_new_mapstd_srvs/EmptyThe node will begin a new map
backupstd_srvs/EmptyBackup the database to "database_path.back" (default ~/.ros/rtabmap.db.back)
set_mode_localizationstd_srvs/EmptySet localization mode
set_mode_mappingstd_srvs/EmptySet mapping mode
set_labelrtabmap_ros/SetLabelSet a label to latest node or a specified node.
set_goalrtabmap_ros/SetGoalSet a topological goal (a node id or a node label in the graph).
octomap_fulloctomap_msgs/GetOctomapGet an OctoMap. Available only if rtabmap_ros is built with octomap.
octomap_binaryoctomap_msgs/GetOctomapGet an OctoMap. Available only if rtabmap_ros is built with octomap.

9.4.4、Parameters

NameTypeDefault valueAnalyze
subscribe_depthbooltrueSubscribe to depth image
subscribe_scanboolfalseSubscribe to laser scan
subscribe_scan_cloudboolfalseSubscribe to laser scan point cloud
subscribe_stereoboolfalseSubscribe to stereo images
subscribe_rgbdboolfalseSubsribe to rgbd_image topic
frame_idstringbase_linkThe frame attached to the mobile base.
map_frame_idstringmapThe frame attached to the map.
odom_frame_idstring‘ ’The frame attached to odometry.
odom_tf_linear_variancedouble0.001When odom_frame_id is used, the first 3 values of the diagonal of the 6x6 covariance matrix are set to this value.
odom_tf_angular_variancedouble0.001When odom_frame_id is used, the last 3 values of the diagonal of the 6x6 covariance matrix are set to this value.
queue_sizeint10Size of message queue for each synchronized topic.
publish_tfbooltruePublish TF from /map to /odom.
tf_delaydouble0.05 
tf_prefixstring‘ ’Prefix to add to generated tf.
wait_for_transformbooltrueWait (maximum wait_for_transform_duration sec) for transform when a tf transform is not still available.
wait_for_transform_durationdouble0.1Wait duration for wait_for_transform.
config_pathstring‘ ’Path of a config files containing RTAB-Map's parameters. Parameters set in the launch file overwrite those in the config file.
database_pathstring.ros/rtabmap.dbPath of the RTAB-Map's database.
gen_scanboolfalseGenerate laser scans from depth images (using the middle horizontal line of the depth image). Not generated if subscribe_scan or subscribe_scan_cloud are true.
gen_scan_max_depthdouble4.0Maximum depth of the laser scans generated.
approx_syncboolfalseUse approximate time synchronization of input messages. If false, note that the odometry input must have also exactly the same timestamps than the input images.
rgbd_camerasint1Number of RGB-D cameras to use (when subscribe_rgbd is true). Well for now, a maximum of 4 cameras can be synchronized at the same time.
use_action_for_goalboolfalseUse actionlib to send the metric goals to move_base.
odom_sensor_syncboolfalseAdjust image and scan poses relatively to odometry pose for each node added to graph.
gen_depthboolfalseGenerate depth image from scan_cloud projection into RGB camera, taking into account displacement of the RGB camera accordingly to odometry and lidar frames.
gen_depth_decimationint1Scale down image size of the camera info received (creating smaller depth image).
gen_depth_fill_holes_sizeint0Fill holes of empty pixels up to this size. Values are interpolated from neighbor depth values. 0 means disabled.
gen_depth_fill_iterationsdouble0.1Maximum depth error (m) to interpolate.
gen_depth_fill_holes_errorint1Number of iterations to fill holes.
map_filter_radiusdouble0.0Filter nodes before creating the maps. Only load data for one node in the filter radius (the latest data is used) up to filter angle (map_filter_angle).
map_filter_angledouble30.0Angle used when filtering nodes before creating the maps. See also map_filter_radius. Used for all published maps.
map_cleanupbooltrueIf there is no subscription to any map cloud_map, grid_map or proj_map, clear the corresponding data.
latchbooltrueIf true, the last message published on the map topics will be saved and sent to new subscribers when they connect.
map_always_updatebooltrueAlways update the occupancy grid map even if the graph has not been updated
map_empty_ray_tracingbooltrueDo ray tracing to fill unknown space for invalid 2D scan's rays (assuming invalid rays to be infinite). Used only when map_always_update is also true.

9.4.5、tf transform

Preparation:

Provide:

map → odom

9.5、Node rtabmapviz

This node starts the visualization interface of RTAB-Map. It is a wrapper for the RTAB-MapGUI library. Its purpose is the same as rviz, but with RTAB-Map specific options.

RGB-D Mapping

9.5.1、Subscribed Topics

NameTypeAnalyze
odomnav_msgs/OdometryOdometry stream. Required if parameters subscribe_depth or subscribe_stereo are true and odom_frame_id is not set.
rgb/imagesensor_msgs/ImageRGB/Mono image. Should be rectified when subscribe_depth is true. Not required if parameter subscribe_stereo is true (use left/image_rect instead).
rgb/camera_infosensor_msgs/CameraInfoRGB camera metadata. Not required if parameter subscribe_stereo is true (use left/camera_info instead).
depth/imagesensor_msgs/ImageRegistered depth image. Required if parameter subscribe_depth is true.
scansensor_msgs/LaserScanLaser scan stream. Required if parameter subscribe_scan is true.
scan_cloudsensor_msgs/PointCloud2Laser scan stream. Required if parameter subscribe_scan_cloud is true.
left/image_rectsensor_msgs/ImageLeft RGB/Mono rectified image. Required if parameter subscribe_stereo is true.
left/camera_infosensor_msgs/CameraInfoLeft camera metadata. Required if parameter subscribe_stereo is true.
right/image_rectsensor_msgs/ImageRight Mono rectified image. Required if parameter subscribe_stereo is true.
right/camera_infosensor_msgs/CameraInfoRight camera metadata. Required if parameter subscribe_stereo is true.
odom_infortabmap_ros/OdomInfoOdometry info. Required if parameter subscribe_odom_info is true.
infortabmap_ros/InfoRTAB-Map's statistics info.
mapDatartabmap_ros/MapDataRTAB-Map's graph and latest node data.
rgbd_imagertabmap_ros/RGBDImageRGB-D synchronized image, only when subscribe_rgbd is true.

9.5.2、Parameters

ParametersTypeDefault valueAnalyze
subscribe_depthboolfalseSubscribe to depth image
subscribe_scanboolfalseSubscribe to laser scan
subscribe_scan_cloudboolfalseSubscribe to laser scan point cloud
subscribe_stereoboolfalseSubscribe to stereo images
subscribe_odom_infoboolfalseSubscribe to odometry info messages
subscribe_rgbdboolfalseSubsribe to rgbd_image topic.
frame_idstringbase_linkThe frame attached to the mobile base.
odom_frame_idstring‘ ’The frame attached to odometry. If empty, rtabmapviz will subscribe to odom topic to get odometry. If set, odometry is got from tf.
tf_prefixstring‘ ’Prefix to add to generated tf.
wait_for_transformboolfalseWait (maximum 1 sec) for transform when a tf transform is not still available.
queue_sizeint10Size of message queue for each synchronized topic.
rgbd_camerasint1Number of RGB-D cameras to use (when subscribe_rgbd is true). Well for now, a maximum of 4 cameras can be synchronized at the same time.

9.5.3、Required tf Transforms